Note: This tutorial assumes that you have completed the previous tutorials: Getting Started with gpsd_client (C++), Beginner Level Tutorials and Publishers and Subscribers. |
Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags. |
Writing a Subscriber for gpsd_client (C++)
Description: This tutorial illustrates a sample code in C++ to get gps data using gpsd_client. We use class methods to bring the gps data to the main function.Tutorial Level: INTERMEDIATE
Contents
Hardware Requirements
This tutorial has been tested with the following devices:
* Garmin 18-18x, 1-5hz LVC (serial connection)
Preliminary Set-Up
Be sure that your GPS is properly connected and working.
Please follow the steps indicated in section 1.5 of Getting Started with gpsd_client (C++).
Creating the Package
Let us start creating a new package for our application called gps_test_pkg which should depend on the package gpsd_client,
$ sudo roscreate-pkg gps_test_pkg gpsd_client
The Code
Now, go to the main folder of the gps_test-pkg package,
$ roscd gps_test_pkg
and create the src folder,
$ mkdir src
Use your favorite text editor to create a file named gpsTest.cpp and copy and paste the following C++ code on it.
// Originally located at: // http://controls.ece.unm.edu/documents/gpsTest.cpp #include <iostream> #include <ros/ros.h> #include <gps_common/GPSFix.h> class GpsTest { public: // Type for GPS messages gps_common::GPSFix gpsMsg; // Constructor GpsTest(ros::NodeHandle nh_) : n(nh_) { // Subscribing to the topic /fix gps_sub = n.subscribe("/fix", 100, &GpsTest::gpsCallback, this); } // Callback Function for the GPS void gpsCallback(const gps_common::GPSFixConstPtr &msg) { gpsMsg = *msg; } private: // Nodehandle ros::NodeHandle n; // Subscriber ros::Subscriber gps_sub; }; int main(int argc, char** argv) { // Variables to store the Latitude and Longitude from the GPS respectively double gpsLat = 0; double gpsLong = 0; // Initializing the node for the GPS ros::init(argc, argv, "gps_Subscriber"); ros::NodeHandle nh_; GpsTest *p = new GpsTest(nh_); // Getting the data from the GPS gpsLong = p->gpsMsg.longitude; gpsLat = p->gpsMsg.latitude; std::cout << "Current Latitude: " << gpsLat << std::endl; std::cout << "Current Longitude " << gpsLong << std::endl; ros::spin(); return 0; }
Compiling the Package
Now, go to the main folder of the package and use your favorite text editor to add the following line to the CMakeList.txt file,
rosbuild_add_executable(gpsTest src/gpsTest.cpp)
Now, proceed to compile the package
$ sudo rosmake --rosdep-install
Running the Node
Now, you should be able to run the node
$ rosrun gps_test_pkg gpsTest
and visualize the latitude and longitude given by the GPS on the terminal.
The Code Explained
Let us put the code in pieces to make it clear.
This section is for including the necessary C++ libraries and packages.
#include <iostream> #include <ros/ros.h> #include <gps_common/GPSFix.h>
In this part of the code we are declaring a class containing all the functions and variables we need to subscribe to the topic containing the GPS data.
class GpsTest {
Here we start declaring the public attributes of the class. The variable gpsMsg stores the GPS data so we can access it from the main function.
public: // Type for GPS messages gps_common::GPSFix gpsMsg;
In this case the constructor of the class is the function which allows us to encapsulate the subscriber gps_sub. We subscribe the node to the /fix topic using a callback of type class method (check section 2.3.2 at Publishers and Subscribers). Since we are encapsulating the node handle n we pass the nodehandle nh_ from the main function via member initializers to the constructor. The colon (:) in the header separates the input parameter from the member initializer.
// Constructor GpsTest(ros::NodeHandle nh_) : n(nh_) { // Subscribing to the topic /fix gps_sub = n.subscribe("/fix", 100, &GpsTest::gpsCallback, this); }
This is the callback signature (check section 2.2 at Publishers and Subscribers) for the callback associated to the GPS. Notice that this callback puts the information data from the GPS in the public variable gpsMsg.
// Callback Function for the GPS void gpsCallback(const gps_common::GPSFixConstPtr &msg) { gpsMsg = *msg; }
We encapsulate the nodehandle n and the subscriber gps_sub by declaring them private variables in the class.
private: // Nodehandle ros::NodeHandle n; // Subscriber ros::Subscriber gps_sub; };
Here is where the main function starts.
int main(int argc, char** argv) {
This section initializes the node with the label gps_Subscriber and declares the nodehandle nh_.
// Initializing the node for the GPS ros::init(argc, argv, "gps_Subscriber"); ros::NodeHandle nh_;
the new operator assigns a storage of the proper size for the object p of type GpsTest by calling the constructor to initialize the object and returning a pointer to the type GpsTest.
GpsTest *p = new GpsTest(nh_);
We use the arrow (->) operator to access the member gpsMsg of the class GpsTest to get the latitude and longitude values from the GPS. We proceed to show the data on the terminal by using the conventional std::cout commands in lines 59 and 60. Finally the ros::spin command waits for new messages from the GPS to run the callback.
// Getting the data from the GPS gpsLong = p->gpsMsg.longitude; gpsLat = p->gpsMsg.latitude; std::cout << "Current Latitude: " << gpsLat << std::endl; std::cout << "Current Longitude " << gpsLong << std::endl; ros::spin(); return 0; }
For a list of the available data given by the gps_common/GPSFix messages besides latitude and longitude, check gps_common/GPSFix.